Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

can: add CAN FD support to STM32G4 and native architecture #20428

Open
wants to merge 9 commits into
base: master
Choose a base branch
from

Conversation

gdoffe
Copy link
Contributor

@gdoffe gdoffe commented Feb 23, 2024

Contribution description

Until now RIOT supports CAN 2.0B. CAN FD increases the payload from 8 to 64 bytes and allows bit rate switching between headers (max. 1Mbits/s) and datas (max. 8Mbits/s).

RIOT supports some architecture featuring CAN FD but there was no drivers for it. That's the case of the STM32G4 family.
Working completely differently than other STM32 featuring CAN 2.0B, I developed a new driver inspired of the existing can driver.

RIOT is aligned on SocketCAN data structures which already handles CAN FD frame, allowing to enable it for native architecture too.

Testing procedure

With nucleo-g431rb board:

# On the nucleo-g431rb
make -C tests/sys/conn_can/ BOARD=nucleo-g431rb -j flash
picocom -b 115200 --imap lfcrlf /dev/ttyACM0

# On a Raspberry Pi4
# Copy attached script test_fdcan.py and follow procedure in comments at the beginning of the script
# Then launch the script
chmod +x test_fdcan.py
./test_fdcan.py

The test_fdcan.py will send a frame with a payload of 64 bytes with the ID 0x77.
On the nucleo-g431rb, start receiving the frame by listening on thread 0, with no timeout:

> test_can recv 0 0 0 77
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F
0: can_stm32_0 77  [40]  00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F

From the nucleo-g431rb, to send a CAN FD frame to the Pi4:

> test_can fdsend 0 10 0 1 2 3 4 5 6 7 8 9 A B C D E F 10 11 12 13 14 15 16 17 18 19 1A 1B 1C 1D 1E 1F 20 21 22 23 24 25 26 27 28 29 2A 2B 2C 2D 2E 2F 30 31 32 33 34 35 36 37 38 39 3A 3B 3C 3D 3E 3F

Output on the Pi4:

$ ./test_fdcan.py 
Python 3.9.2
Press CTL-C to exit

Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]
 Rx 0x40 bytes with ID=0x10 is_fd=True: 0x0 0x1 0x2 0x3 0x4 0x5 0x6 0x7 0x8 0x9 0xa 0xb 0xc 0xd 0xe 0xf 0x10 0x11 0x12 0x13 0x14 0x15 0x16 0x17 0x18 0x19 0x1a 0x1b 0x1c 0x1d 0x1e 0x1f 0x20 0x21 0x22 0x23 0x24 0x25 0x26 0x27 0x28 0x29 0x2a 0x2b 0x2c 0x2d 0x2e 0x2f 0x30 0x31 0x32 0x33 0x34 0x35 0x36 0x37 0x38 0x39 0x3a 0x3b 0x3c 0x3d 0x3e 0x3f 
Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]
Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]
Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]
Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]
Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]
Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]
Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]
Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]
 Rx 0x40 bytes with ID=0x10 is_fd=True: 0x0 0x1 0x2 0x3 0x4 0x5 0x6 0x7 0x8 0x9 0xa 0xb 0xc 0xd 0xe 0xf 0x10 0x11 0x12 0x13 0x14 0x15 0x16 0x17 0x18 0x19 0x1a 0x1b 0x1c 0x1d 0x1e 0x1f 0x20 0x21 0x22 0x23 0x24 0x25 0x26 0x27 0x28 0x29 0x2a 0x2b 0x2c 0x2d 0x2e 0x2f 0x30 0x31 0x32 0x33 0x34 0x35 0x36 0x37 0x38 0x39 0x3a 0x3b 0x3c 0x3d 0x3e 0x3f 
Message sent ID=0x77, Datas=[0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63]

On the native architecture, you can reproduce the same test by setting up virtual can interface:

#!/bin/bash                                                                     
                                                                                
# vcan0                                                                         
sudo ip link delete vcan0                                                       
# To bring up CAN FD interface mtu size must increased to 72                    
sudo ip link add dev vcan0 type vcan bitrate 500000 dbitrate 1000000 fd on sample-point 0.875 mtu 72 
sudo ip link set up vcan0 

test_fdcan.py.zip

@github-actions github-actions bot added Platform: native Platform: This PR/issue effects the native platform Platform: ARM Platform: This PR/issue effects ARM-based platforms Area: tests Area: tests and testing framework Area: build system Area: Build system Area: drivers Area: Device drivers Area: boards Area: Board ports Platform: ESP Platform: This PR/issue effects ESP-based platforms Area: cpu Area: CPU/MCU ports Area: sys Area: System Area: Kconfig Area: Kconfig integration labels Feb 23, 2024
@gdoffe gdoffe changed the title Add CAN FD support to STM32G4 and native architecture can: add CAN FD support to STM32G4 and native architecture Feb 23, 2024
@benpicco benpicco requested a review from wosym February 27, 2024 09:58
canid_t can_id; /**< 32 bit CAN_ID + EFF/RTR/ERR flags */
uint8_t can_dlc; /**< frame payload length in byte (0 .. CAN_MAX_DLEN) */
uint8_t len; /**< frame payload length in byte (0 .. CAN_MAX_DLEN) */
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why not keep it dlc and have a function that calculate len from dlc and backward

this change requires all users and drivers to change

Copy link
Contributor

@kfessel kfessel Mar 8, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

https://www.kernel.org/doc/html/latest/networking/can.html

seems like they went with a union and a separate fd_canframe type

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Because as I explain in my commit message, can_dlc is deprecated. It is explained also inside the link you provide:

Remark: The len element contains the payload length in bytes and should be used instead of can_dlc.
The deprecated can_dlc was misleadingly named as it always contained the plain payload length
in bytes and not the so called 'data length code' (DLC).

My first commit already does that change from can_dlc to len for whole RIOT components.
It then allows native architecture to use canfd_frame from libsocketcan which does not allow deprecated can_dlc.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

'struct can_frame' is not deprecated ( and it still contains the dlc field ( that one is deprecated) (in union to len))
socket can has a new separate struct canfd_frame that does not replace struct can_frame.

esspecially on embedded systems its a good idea to keep separate lean structure definitions around. (every canfd_fame you prepare takes 64 + 8 bytes while a can_frame only takes 16 if you need some can_fd messages but many can_messages there will be a huge amount of "wasted" memory"

there are messages that one just might want to keep around and not generate:
switch motor on 16 bytes or 72 bytes
switch motor off 16 bytes or 72 bytes
emegency stop 16 bytes or 72 bytes
...

before this PR on can have a "struct can_frame" that is working on linux and use it on RIOT

after this pr "struct can_frame" is not available if "MODULE_FDCAN" is active

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good catch, I fixed the PR in this way, being able to use struct can_frame when fdcan module is enabled.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

now the user can access struct can_frame but they wont be able to use it because every function is still expecting struct canfd_frame ( through the typedef)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As SocketCAN documentaion (till the link you mentioned before) says:

The struct canfd_frame and the existing struct can_frame have the can_id, the payload length and the
payload data at the same offset inside their structures. This allows to handle the different
structures very similar. When the content of a struct can_frame is copied into a struct canfd_frame
all structure elements can be used as-is - only the data[] becomes extended.

So a user can use a struct can_frame at the price of a cast to can_frame_t or struct canfd_frame.

The documentation also says:

When introducing the struct canfd_frame it turned out that the data length code (DLC) of the
struct can_frame was used as a length information as the length and the DLC has a 1:1 mapping
in the range of 0 .. 8. To preserve the easy handling of the length information the canfd_frame.len
element contains a plain length value from 0 .. 64. So both canfd_frame.len and can_frame.len
are equal and contain a length information and no DLC.

So the only risk would be to have a len upper than 8 for a struct can_frame but the risk is reasonable as it should be handled by the driver. It was not the case for this PR but just added a fixup commit for this 😅

(I will test it in couple of days as I do not have my nucleo-g431rb now).

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So i was able to test sending struct can_frame by modifying tests/sys/conn_can/main.c in that way:

diff --git a/tests/sys/conn_can/main.c b/tests/sys/conn_can/main.c
index b470a63689..3712c697dc 100644
--- a/tests/sys/conn_can/main.c
+++ b/tests/sys/conn_can/main.c
@@ -138,7 +138,8 @@ static int _send(int argc, char **argv, bool rtr)
         print_usage();
         return 1;
     }
-    can_frame_t frame;
+    struct can_frame frame = { 0 };
+
     int ifnum = strtol(argv[2], NULL, 0);
     if (ifnum >= CAN_DLL_NUMOF) {
         puts("Invalid interface number");
@@ -152,7 +153,7 @@ static int _send(int argc, char **argv, bool rtr)
         frame.can_id = strtoul(argv[3], NULL, 16);
         frame.len = argc - 4;
     }
-    if (frame.len > DEFAULT_CAN_MAX_DLEN) {
+    if (frame.len > CAN_MAX_DLEN) {
         puts("Invalid length");
         return 1;
     }
@@ -166,13 +167,10 @@ static int _send(int argc, char **argv, bool rtr)
             frame.data[i] = strtol(argv[4 + i], NULL, 16);
         }
     }
-#ifdef MODULE_FDCAN
-    frame.flags |= CANFD_BRS | CANFD_FDF;
-#endif
 
     conn_can_raw_t conn;
     conn_can_raw_create(&conn, NULL, 0, ifnum, 0);
-    int ret = conn_can_raw_send(&conn, &frame, 0);
+    int ret = conn_can_raw_send(&conn, (can_frame_t*)&frame, 0);
     if (ret < 0) {
         puts("Error when trying to send");
     }

On the nucleo:

> test_can send 0 10 20 30

On the Pi4:

Rx 0x2 bytes with ID=0x10 is_fd=False: 0x20 0x30

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

My first commit already does that change from can_dlc to len for whole RIOT components.
It then allows native architecture to use canfd_frame from libsocketcan which does not allow deprecated can_dlc.

  • but it doesn't do that in users application
  • it does not change hunderts of books written about classic can its frames
  • code that just needs classic can
    and there dlc is the name for the field that contains the number of bytes (up to 8).

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done

Comment on lines 731 to 742
can->NBTP &= ~FDCAN_NBTP_NSJW;
can->NBTP |= (dev->candev.bittiming.sjw - 1) << FDCAN_NBTP_NSJW_Pos;
/* Phase Seg 2 */
can->NBTP &= ~FDCAN_NBTP_NTSEG2;
can->NBTP |= (dev->candev.bittiming.phase_seg2 - 1) << FDCAN_NBTP_NTSEG2_Pos;
/* Phase Seg 1 */
can->NBTP &= ~FDCAN_NBTP_NTSEG1;
can->NBTP |= (dev->candev.bittiming.phase_seg1
+ dev->candev.bittiming.prop_seg - 1) << FDCAN_NBTP_NTSEG1_Pos;
/* BRP */
can->NBTP &= ~FDCAN_NBTP_NBRP;
can->NBTP |= (dev->candev.bittiming.brp - 1) << FDCAN_NBTP_NBRP_Pos;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

multiple writes can be avoided here

and for the other registers as well

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done

__func__, get_channel_id(can), can->TDCR);
}

static uint32_t fddlc_to_dlc(__uint32_t fddlc) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

if dlc is wrong in the struct can_frame it is even more wrong in this function name, i mean it is not dlc that is wrong but fddlc since that is len while dlc is dlc the dlc of a fd frame does not represent its len

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

static functions in riot usually strat with an _

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

if dlc is wrong in the struct can_frame it is even more wrong in this function name, i mean it is not dlc that is wrong but fddlc since that is len while dlc is dlc the dlc of a fd frame does not represent its len

Completly right, I noticed that after the last push, already fixed it but not pushed yet, I will do it with other fixes.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done

@kfessel kfessel added the Process: API change Integration Process: PR contains or issue proposes an API change. Should be handled with care. label Mar 21, 2024
@gdoffe gdoffe requested a review from kfessel March 23, 2024 00:30
frame.data[i] = strtol(argv[4 + i], NULL, 16);
}
}
#ifdef MODULE_FDCAN
frame.flags |= CANFD_BRS | CANFD_FDF;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this test should be able to send non FD frames even if the hardware supports fd frames

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

on a short look 44.3.2 of the manual seems to me like enabling these bits will transfer the frame in fd mode -> this function only sends fd frames if the module_fdcan is used

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That's correct, thus that means that if you want to send non FD frames when MODULE_FDCAN is used, you cannot (as you mention in your previous answer).

My first idea is to add an option to command test_can send to choose between for FD or non FD frame.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe add a new function that sends fd frames and let the old one send can-classic frames

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

eg test_can send test_can fdsend they can both be hadled by the send function which decides by string matching whether to set or not set the fd flags

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ok, seems good to me.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done.:)

@benpicco benpicco added the CI: ready for build If set, CI server will compile all applications for all available boards for the labeled PR label Mar 27, 2024
@riot-ci
Copy link

riot-ci commented Mar 27, 2024

Murdock results

✔️ PASSED

3347170 tests/conn_can: make test support CAN FD

Success Failures Total Runtime
10215 0 10215 19m:21s

Artifacts

@gdoffe
Copy link
Contributor Author

gdoffe commented Apr 9, 2024

I noticed some problems around filtering, not sure where it comes from, I have to check. But just to inform it is not full ready yet.

@benpicco
Copy link
Contributor

I noticed some problems around filtering, not sure where it comes from, I have to check.

Any news on that? 🙂

@gdoffe
Copy link
Contributor Author

gdoffe commented Oct 8, 2024

I noticed some problems around filtering, not sure where it comes from, I have to check.

Any news on that? 🙂

Yes. Filters management got bugs, I had to rewrite it.

main problem was the management of standard and extended filters and also the default policy when no filters applied to the incoming frames. Non matching frames were accepted, instead of rejected.

It is fixed now.

I also modified the test to automatically add an "accept all frames" filter when no filters is specified:
image

In this screenshot, as you can see, first thread is receiving all CAN frames and second thread only those with ID 0x10000.

Displaying filters is working also:

> test_can get_filter 0
Filter 0: 0x0
Mask 0: 0x0
Filter 1: 0x10000
Mask 1: 0x1fffffff

When I close the receiving thread, filters are well removed:

> test_can close 0
0: recv terminated: ret=-113
> test_can get_filter 0
Filter 0: 0x10000
Mask 0: 0x1fffffff

"Reactivating" the receiving thread creates a filter again:

> test_can recv 0 0 0 77 78 79 80
> test_can get_filter 0
Filter 0: 0x77
Mask 0: 0x7ff
Filter 1: 0x78
Mask 1: 0x7ff
Filter 2: 0x79
Mask 2: 0x7ff
Filter 3: 0x80
Mask 3: 0x7ff
Filter 4: 0x10000
Mask 4: 0x1fffffff

Closing the receiving thread again deletes all its related filters:

> test_can close 0
0: recv terminated: ret=-113
> test_can get_filter 0
Filter 0: 0x10000
Mask 0: 0x1fffffff

@gdoffe
Copy link
Contributor Author

gdoffe commented Oct 8, 2024

An other concern is the mandatory hardware parameter that cannot have a default value CONFIG_FDCAN_DEVICE_TRANSCEIVER_LOOP_DELAY.

I force it to a fake value of 0 when in CI to avoid undefined macro when tests build (when RIOT_CI_BUILD is set to 1).

However, I did the setup of this variable through Kconfig also and I do not know if it the best way to do it.

@gdoffe gdoffe requested a review from kfessel October 22, 2024 21:42
gdoffe and others added 9 commits November 3, 2024 22:16
RIOT implementation of CAN bus relies on SocketCAN model.
Since commit c398e56 (can: add optional DLC element to Classical CAN
frame structure), '__u8 can_dlc' attribute of struct can_frame is
considered as deprecated in SocketCAN and kept for legacy support.
Attribute '__u8 len' should be used instead.

	union {
		/* CAN frame payload length in byte (0 .. CAN_MAX_DLEN)
		 * was previously named can_dlc so we need to carry that
		 * name for legacy support
		 */
		__u8 len;
		__u8 can_dlc; /* deprecated */
	};

Moreover, CAN FD frame structure does not support legacy attribute
'can_dlc', making 'len' mandatory for incoming CAN FD support in RIOT.

	struct canfd_frame {
		canid_t can_id;  /* 32 bit CAN_ID + EFF/RTR/ERR flags */
		__u8    len;     /* frame payload length in byte */
		__u8    flags;   /* additional flags for CAN FD */
		__u8    __res0;  /* reserved / padding */
		__u8    __res1;  /* reserved / padding */
		__u8    data[CANFD_MAX_DLEN]
__attribute__((aligned(8)));
	};

Signed-off-by: Gilles DOFFE <[email protected]>
Whole CAN code in RIOT is using 'struct can_frame' to represent a CAN
frame.
However incoming CAN FD support will bring 'struct canfd_frame' to
represent CAN FD frames.
Even if the 'struct canfd_frame' has additional flags and a bigger
payload, it is aligned on 'struct can_frame' and thus they can be
referenced by the same pointers in the code.

As it is impossible to predict which one will be used in RIOT, just
define a new type 'can_frame_t' which will map to the right struct
according to the MCU CAN supported format.

Signed-off-by: Gilles DOFFE <[email protected]>
This pseudomodule is used to enable code depending on CAN FD support.

Signed-off-by: Gilles DOFFE <[email protected]>
Add CAN FD specifities to CAN system library in RIOT:
* 64 bytes payload
* Bit rate switching
* Error State Indicator

Signed-off-by: Gilles DOFFE <[email protected]>
During the data phase of a FDCAN transmission only one node is
transmitting, all others are receivers. The length of the bus line has
no impact.
When transmitting via pin FDCAN_TX the protocol controller receives the
transmitted data from its local CAN transceiver via pin FDCAN_RX. The
received data is delayed by the CAN transceiver loop delay.
If this delay is greater than TSEG1 (time segment before sample point),
a bit error is detected. Without transceiver delay compensation, the bit
rate in the data phase of a FDCAN frame is limited by the transceiver's
loop delay.

Since this parameter is related to the transceiver used, there cannot be
a default value, and it must be explicitly defined with the
configuration variable CONFIG_FDCAN_DEVICE_TRANSCEIVER_LOOP_DELAY.

Signed-off-by: Gilles DOFFE <[email protected]>
Until now, STM32 MCUs classic CAN support is coded in can.c file.
However CAN FD in STM32G4 family is designed in a very different way:
* CAN FD channels are independant
* CAN FD channel configuration is done in a dedicated RAM block called
  message RAM, with one message RAM per channel
* Each message RAM is divided this way:
  - 11-bit filter (28 elements / 28 words)
  - 29-bit filter (8 elements / 16 words)
  - Rx FIFO 0 (3 elements / 54 words)
  - Rx FIFO 1 (3 elements / 54 words)
  - Tx event FIFO (3 elements / 6 words)
  - Tx buffers (3 elements / 54 words)

Due to these design differences with other STM32 MCUs, the choice is
made to split the driver in two files:
* classiccan.c for STM32 MCUs that support classical CAN. This file
  has just been renamed (previously can.c) to avoid build conflicts
  but does not introduce changes
* fdcan.c for STM32 MCUs that support CAN FD

Message RAM definitions is not provided in CMSIS headers of the STM32G4
family, they are defined in fdcandev_stm32.h. Those definitions could be
extracted to a new file for each STM32 families as some differences
exist with other STM32 families that support CAN FD (for instance
STM32H7). This could be done in a futher commit, according to new
families requirements.

CAN hardware parameters stay similar and are kept in can_params.h.

There are 36 filters per channel:
* 28 first filters are standard ID (11 bit) filters
* 8 last filters are extended ID (29 bit) filters

On each Tx frame sent, the STM32G4 can store Tx events in a dedicated
FIFO. This feature is not yet implemented and Tx event FIFO is disabled
by default.
Automatic retransmission on arbitration loss is enabled by default by
the STM32G4.

About Rx, if no filter is configured, all frames are accepted by
default.

Signed-off-by: Gilles DOFFE <[email protected]>
As CAN FD is already supported by SocketCAN on Linux, just enable the
fdcan pseudomodule and allow CAN FD frames.

Signed-off-by: Gilles DOFFE <[email protected]>
Enable periph_can to add CAN FD support to nucleo-g431rb.

Signed-off-by: Gilles DOFFE <[email protected]>
Increase Shell buffer size for 64 bytes payload length of CAN FD frame.
This also implies to increase main thread stack size and especially for
native architectures.
Add two new sub-commands to test_can command:
* fdsend: to send a CAN FD frame
* fdsendrtr: to send a CAN FD RTR frame (payload length = 0).

Signed-off-by: Gilles DOFFE <[email protected]>
@gdoffe
Copy link
Contributor Author

gdoffe commented Nov 5, 2024

I squashed every thing here, so on my side thats ready to be merged. 😉

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Area: boards Area: Board ports Area: build system Area: Build system Area: cpu Area: CPU/MCU ports Area: drivers Area: Device drivers Area: Kconfig Area: Kconfig integration Area: sys Area: System Area: tests Area: tests and testing framework CI: ready for build If set, CI server will compile all applications for all available boards for the labeled PR Platform: ARM Platform: This PR/issue effects ARM-based platforms Platform: ESP Platform: This PR/issue effects ESP-based platforms Platform: native Platform: This PR/issue effects the native platform Process: API change Integration Process: PR contains or issue proposes an API change. Should be handled with care.
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants